In [1]:
using AutomotiveDrivingModels
using AutoViz
using EzXML
using AutoUrban
WARNING: Method definition copy!(Array{Float64, 1}, AutomotiveDrivingModels.LatLonAccel) in module AutomotiveDrivingModels at /home/eric/.julia/v0.6/AutomotiveDrivingModels/src/2d/actions/lat_lon_accel.jl:13 overwritten in module AutoUrban at /home/eric/.julia/v0.6/AutoUrban/src/simulation/actions.jl:10.
In [2]:
#Add segments
roadway = Roadway()
origin = VecSE2(-50.0,0.0,0.0)
laneLength = 30.0
nlanes = 4
add_line!(origin,nlanes,laneLength,roadway)
origin = VecSE2(0.0,-20.0,-0.4*pi)
laneLength = 30.0
nlanes = 4
add_line!(origin,nlanes,laneLength,roadway)
origin = VecSE2(15.0,8.0,0.2*pi)
laneLength = 30.0
nlanes = 4
add_line!(origin,nlanes,laneLength,roadway)
origin = VecSE2(5.0,20.0,0.4*pi)
laneLength = 30.0
nlanes = 4
add_line!(origin,nlanes,laneLength,roadway)
roadway
Out[2]:
In [3]:
#Specify connections
#A Junction contains several Connections
#Connection(1,3) means connect all lanes from segment 1 to segment 3
#Connection(1,2,0,[(1,1),(2,2)]) means connect segment 1 and 2 from lane 1 in segment 1 to lane 2 in segment 2,
#lane 2 in segment 1 to lane 2 in segment2
junctions=[Junction([Connection(1,2,0,[(1,1),(2,2)]),Connection(1,3),Connection(1,4)])]
Out[3]:
1-element Array{AutoUrban.Junction,1}:
AutoUrban.Junction(AutoUrban.Connection[AutoUrban.Connection(1, 2, 0, Tuple{Int64,Int64}[(1, 1), (2, 2)]), AutoUrban.Connection(1, 3, 0, Tuple{Int64,Int64}[]), AutoUrban.Connection(1, 4, 0, Tuple{Int64,Int64}[])])
In [4]:
#Add all junctions
for junction in junctions
add_junction!(junction,roadway)
end
roadway
Out[4]:
In [5]:
#Initialze
doc,r = initialize_XML()
#Convert roadway and ignoring any junctions
convert_roadway!(r,roadway)
#Handle junctions
handle_junctions(r,junctions,roadway)
prettyprint(doc)
<?xml version="1.0" encoding="UTF-8"?>
<OpenDRIVE>
<header revMajor="1" revMinor="4" name="" version="1.00" data="Tue Mar 21 15:00:43 2017" north="0" south="0" east="0" west="0"></header>
<road name="" id="1" length="30.0" junction="-1">
<type s="0" type="rural"/>
<link><successor elementType="junction" elementId="1"/></link>
<planView>
<geometry s="0.0" x="-50.0" y="0.0" hdg="0.0" length="30.0">
<line/>
</geometry>
</planView>
<lanes>
<laneOffset s="0.0" a="10.5" b="0" c="0" d="0"/>
<laneSection s="0">
<left/>
<center>
<lane id="0" type="driving" level="false"><roadMark sOffset="0.0" type="solid" weight="standard" color="standard" width="0.5" laneChange="both"/></lane>
</center>
<right>
<lane id="-4" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link></link>
</lane>
<lane id="-3" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link></link>
</lane>
<lane id="-2" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link></link>
</lane>
<lane id="-1" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link></link>
</lane>
</right>
</laneSection>
</lanes>
</road>
<road name="" id="2" length="30.0" junction="-1">
<type s="0" type="rural"/>
<link><predecessor elementType="road" elementId="6" contactPoint="end"/></link>
<planView>
<geometry s="0.0" x="0.0" y="-20.0" hdg="5.026548245743669" length="30.0">
<line/>
</geometry>
</planView>
<lanes>
<laneOffset s="0.0" a="10.5" b="0" c="0" d="0"/>
<laneSection s="0">
<left/>
<center>
<lane id="0" type="driving" level="false"><roadMark sOffset="0.0" type="solid" weight="standard" color="standard" width="0.5" laneChange="both"/></lane>
</center>
<right>
<lane id="-4" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-2"/></link>
</lane>
<lane id="-3" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-1"/></link>
</lane>
<lane id="-2" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link></link>
</lane>
<lane id="-1" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link></link>
</lane>
</right>
</laneSection>
</lanes>
</road>
<road name="" id="3" length="30.0" junction="-1">
<type s="0" type="rural"/>
<link><predecessor elementType="road" elementId="8" contactPoint="end"/></link>
<planView>
<geometry s="0.0" x="15.0" y="8.0" hdg="0.6283185307179586" length="30.0">
<line/>
</geometry>
</planView>
<lanes>
<laneOffset s="0.0" a="10.5" b="0" c="0" d="0"/>
<laneSection s="0">
<left/>
<center>
<lane id="0" type="driving" level="false"><roadMark sOffset="0.0" type="solid" weight="standard" color="standard" width="0.5" laneChange="both"/></lane>
</center>
<right>
<lane id="-4" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-4"/></link>
</lane>
<lane id="-3" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-3"/></link>
</lane>
<lane id="-2" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-2"/></link>
</lane>
<lane id="-1" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-1"/></link>
</lane>
</right>
</laneSection>
</lanes>
</road>
<road name="" id="4" length="30.0" junction="-1">
<type s="0" type="rural"/>
<link><predecessor elementType="road" elementId="10" contactPoint="end"/></link>
<planView>
<geometry s="0.0" x="5.0" y="20.0" hdg="1.2566370614359172" length="30.0">
<line/>
</geometry>
</planView>
<lanes>
<laneOffset s="0.0" a="10.5" b="0" c="0" d="0"/>
<laneSection s="0">
<left/>
<center>
<lane id="0" type="driving" level="false"><roadMark sOffset="0.0" type="solid" weight="standard" color="standard" width="0.5" laneChange="both"/></lane>
</center>
<right>
<lane id="-4" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-4"/></link>
</lane>
<lane id="-3" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-3"/></link>
</lane>
<lane id="-2" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-2"/></link>
</lane>
<lane id="-1" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-1"/></link>
</lane>
</right>
</laneSection>
</lanes>
</road>
<road name="" id="5" length="23.35254706942323" junction="1">
<type s="0" type="rural"/>
<link><predecessor elementType="road" elementId="1" contactPoint="end"/><successor elementType="road" elementId="6" contactPoint="start"/></link>
<planView>
<geometry s="0.0" x="-20.0" y="-3.552713678800501e-15" hdg="0.0" length="23.35254706942323">
<arc curvature="-0.05381156315412381"/>
</geometry>
</planView>
<lanes>
<laneOffset s="0.0" a="4.5" b="0" c="0" d="0"/>
<laneSection s="0">
<left/>
<center>
<lane id="0" type="driving" level="false"><roadMark sOffset="0.0" type="solid" weight="standard" color="standard" width="0.5" laneChange="both"/></lane>
</center>
<right>
<lane id="-2" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-4"/><successor id="-1"/></link>
</lane>
<lane id="-1" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-3"/><successor id="-1"/></link>
</lane>
</right>
</laneSection>
</lanes>
</road>
<road name="" id="6" length="7.527638409423471" junction="-1">
<type s="0" type="rural"/>
<link><predecessor elementType="junction" elementId="1"/><successor elementType="road" elementId="2" contactPoint="start"/></link>
<planView>
<geometry s="0.0" x="-2.326168196021451" y="-12.840790438404124" hdg="5.026548245743669" length="7.527638409423471">
<line/>
</geometry>
</planView>
<lanes>
<laneOffset s="0.0" a="4.5" b="0" c="0" d="0"/>
<laneSection s="0">
<left/>
<center>
<lane id="0" type="driving" level="false"><roadMark sOffset="0.0" type="solid" weight="standard" color="standard" width="0.5" laneChange="both"/></lane>
</center>
<right>
<lane id="-2" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><successor id="-4"/></link>
</lane>
<lane id="-1" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><successor id="-3"/></link>
</lane>
</right>
</laneSection>
</lanes>
</road>
<road name="" id="7" length="10.37853170259797" junction="1">
<type s="0" type="rural"/>
<link><predecessor elementType="road" elementId="1" contactPoint="end"/><successor elementType="road" elementId="8" contactPoint="start"/></link>
<planView>
<geometry s="0.0" x="-20.0" y="0.0" hdg="0.0" length="10.37853170259797">
<line/>
</geometry>
</planView>
<lanes>
<laneOffset s="0.0" a="10.5" b="0" c="0" d="0"/>
<laneSection s="0">
<left/>
<center>
<lane id="0" type="driving" level="false"><roadMark sOffset="0.0" type="solid" weight="standard" color="standard" width="0.5" laneChange="both"/></lane>
</center>
<right>
<lane id="-4" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-4"/><successor id="-1"/></link>
</lane>
<lane id="-3" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-3"/><successor id="-3"/></link>
</lane>
<lane id="-2" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-2"/><successor id="-2"/></link>
</lane>
<lane id="-1" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-1"/><successor id="-1"/></link>
</lane>
</right>
</laneSection>
</lanes>
</road>
<road name="" id="8" length="26.319348306896174" junction="-1">
<type s="0" type="rural"/>
<link><predecessor elementType="junction" elementId="1"/><successor elementType="road" elementId="3" contactPoint="start"/></link>
<planView>
<geometry s="0.0" x="-9.621468297402028" y="0.0" hdg="0.0" length="26.319348306896174">
<arc curvature="0.02387287570313157"/>
</geometry>
</planView>
<lanes>
<laneOffset s="0.0" a="10.5" b="0" c="0" d="0"/>
<laneSection s="0">
<left/>
<center>
<lane id="0" type="driving" level="false"><roadMark sOffset="0.0" type="solid" weight="standard" color="standard" width="0.5" laneChange="both"/></lane>
</center>
<right>
<lane id="-4" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><successor id="-4"/></link>
</lane>
<lane id="-3" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><successor id="-3"/></link>
</lane>
<lane id="-2" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><successor id="-2"/></link>
</lane>
<lane id="-1" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><successor id="-1"/></link>
</lane>
</right>
</laneSection>
</lanes>
</road>
<road name="" id="9" length="32.00060972919534" junction="1">
<type s="0" type="rural"/>
<link><predecessor elementType="road" elementId="1" contactPoint="end"/><successor elementType="road" elementId="10" contactPoint="start"/></link>
<planView>
<geometry s="0.0" x="-20.0" y="0.0" hdg="0.0" length="32.00060972919534">
<arc curvature="0.03926915993383216"/>
</geometry>
</planView>
<lanes>
<laneOffset s="0.0" a="10.5" b="0" c="0" d="0"/>
<laneSection s="0">
<left/>
<center>
<lane id="0" type="driving" level="false"><roadMark sOffset="0.0" type="solid" weight="standard" color="standard" width="0.5" laneChange="both"/></lane>
</center>
<right>
<lane id="-4" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-4"/><successor id="-1"/></link>
</lane>
<lane id="-3" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-3"/><successor id="-3"/></link>
</lane>
<lane id="-2" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-2"/><successor id="-2"/></link>
</lane>
<lane id="-1" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><predecessor id="-1"/><successor id="-1"/></link>
</lane>
</right>
</laneSection>
</lanes>
</road>
<road name="" id="10" length="2.5276384094234707" junction="-1">
<type s="0" type="rural"/>
<link><predecessor elementType="junction" elementId="1"/><successor elementType="road" elementId="4" contactPoint="start"/></link>
<planView>
<geometry s="0.0" x="4.218916775853286" y="17.596073019879892" hdg="1.2566370614359172" length="2.5276384094234707">
<line/>
</geometry>
</planView>
<lanes>
<laneOffset s="0.0" a="10.5" b="0" c="0" d="0"/>
<laneSection s="0">
<left/>
<center>
<lane id="0" type="driving" level="false"><roadMark sOffset="0.0" type="solid" weight="standard" color="standard" width="0.5" laneChange="both"/></lane>
</center>
<right>
<lane id="-4" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><successor id="-4"/></link>
</lane>
<lane id="-3" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><successor id="-3"/></link>
</lane>
<lane id="-2" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><successor id="-2"/></link>
</lane>
<lane id="-1" type="driving" level="false">
<width sOffset="0" a="3.0" b="0.0" c="0.0" d="0.0"/>
<roadMark sOffset="0.0" type="broken" weight="standard" color="standard" width="0.5" laneChange="both"/>
<link><successor id="-1"/></link>
</lane>
</right>
</laneSection>
</lanes>
</road>
<junction name="" id="1">
<connection id="0" incomingRoad="1" connectingRoad="5" contactPoint="start">
<laneLink from="-4" to="-2"/>
<laneLink from="-3" to="-1"/>
</connection>
<connection id="1" incomingRoad="1" connectingRoad="7" contactPoint="start">
<laneLink from="-4" to="-4"/>
<laneLink from="-3" to="-3"/>
<laneLink from="-2" to="-2"/>
<laneLink from="-1" to="-1"/>
</connection>
<connection id="2" incomingRoad="1" connectingRoad="9" contactPoint="start">
<laneLink from="-4" to="-4"/>
<laneLink from="-3" to="-3"/>
<laneLink from="-2" to="-2"/>
<laneLink from="-1" to="-1"/>
</connection>
</junction>
</OpenDRIVE>
In [6]:
#Write out the file
write("test_out.xodr",doc)
Out[6]:
15731
In [ ]:
Content source: sisl/VirtualTestDrive.jl
Similar notebooks: